Skip to content


tag  jupyter  tips  ai  deep learning  beginner  regression  reinforcement learning  q learning  gym  gymnasium  ardupilot  None  ros2  dds  micro ros  xrce  sitl  plugin  SITL  debug  rangefinder  pymavlink  mavros  gazebo  distance sensor  system_time  timesync  cmake  gtest  ctest  101  cpp  c++  format  fmt  multithreading  spdlog  cyclonedds  eprosima  fastdds  simulation  config  ignition  bridge  sdf  ign-transport  camera  sensors  lidar  aptly  apt  repository  repo  local  mirror  encryption  pgp  docker  container  state  networking  network  nvidia  python  app  devcontainer  gui  tutorial  volume  mount  compose  multi-stage  stage  docker compose  git  bundle  submodules  github  hooks  pre-commit  lxd  lxc  x11  profile  vscode  marpit  presentation  marp  markdown  mermaid  mkdocs  video  ffmpeg  gstreamer  cheat-sheet  sdp  v4l2loopback  gi  kml  geo  gis  spatial  gdal  ogr  raster  vector  snippets  cheat Sheet  asyncio  future  click  cli  dev container  deb  debian  package  setup  stdeb  project  hydra  yaml  configuration  numpy  template  black  isort  templates  cookiecutter  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  from a-z  logging  pytest.ini  mock  enum  flag  iterator  generator  yml  logging config  tuple  namedtuple  typing  annotation  generic  literal  protocol  self  typed dict  typevar  pyzmq  zmq  msgpack  action  namespace  remap  control2  ros2_control  effort  velocity  gdb  qos  plugins  msg  node  zero-copy  shm  algorithm  calibration  diff  pid  dev  colcon  colcon_cd  settings  behavior  py_trees  bt  behavior_trees  blackboard  plot  visualization  debugging  diagnostic  DiagnosticTask  diagnostics  tutorials  gst  math  apm  rat_runtime_monitor  bag  rosbag  rosbags  tools  ros  web  rosbridge  vue  binding  discovery  gazebo-classic  launch  spawn  model  cook  gps  imu  ray  gazebo_ros_ray_sensor  ultrsonic  range  ultrasonic  gazebo classic  wrench  odom  ign  gz  xacro  ros_ign  diff_drive  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  nav  slam  test  rclpy  goal abort  cancel goal  action client  action server  custom messages  executor  MultiThreadedExecutor  SingleThreadedExecutor  param  dynamic-reconfigure  service  client  setup.py  package.xml  parameter  parameters  custom  msgs  executers  pub  sub  rqt  rviz  rviz2  pose  marker  tf2  local_setup  rosdep  package manager  project settings  vcstool  urdf  robot_state_publisher  urdf_to_graphiz  joint  link  zenoh  tags  hands on  webinar  cross-compiler  nano  rpi  texture  joints  tmuxp  loop device  rootfs  embedded  zah  linux  rm  ubuntu  sudo  sudoers  nopasswd  visudo  udev  key  gpg  sign  commands  update-alternative  dpkg  ip  ss  netstat  snap  deploy  ssh  systemd  socat  serial  udp  tc  mtu  select  robotics  path planning  trajectory  speed  kalman_filter  kalman  filter  control  code  extensions  json  schema  yocto  poky  qemu  projects  courses to follow  drone  quad  uav  design  vrx  buoyancy 

Part8 - QoS

ROS2 QoS allows users to fine-tune the transmission behavior according to their own applications


Topics in ROS2 have three dimensions:

  • Name: string
  • Type: msg type like std_msgs/String
  • QoS: Define extra promises about the pub/sub behavior

QoS#

  • QoS Policy: QoS “type” or “setting”
  • QoS Profile: A complete group of all policies
  • QoS Offer:
  • QoS Request:
  • Compatibility:
check topic qos settings
ros2 topic info --verbose </topic name>

Policy#

Policy Description
History Keep last: only store up to N samples, configurable via the queue depth option.
Keep all: store all samples, subject to the configured resource limits of the underlying middleware.
Depth Depth of history queue when specifying Keep last
Reliability Best effort: attempt to deliver samples, but may lose them if the network is not robust.
Reliable: guarantee that samples are delivered, may retry multiple times.
Durability Transient local: the publisher becomes responsible for persisting samples for “late-joining” subscribers.
Volatile: no attempt is made to persist samples.
Deadline Duration: the expected maximum amount of time between subsequent messages being published to a topic
Lifespan how long the sent message can live
Liveliness Liveliness sets the Lease Duration, and the publisher is considered offline after a certain time
Automatic
Manual by topic

Profile#

A QoS profile defines a set of policies that are expected to go well together for a particular use case.
for example:

  • service_default
  • sensor_data
  • parameters
  • system_default

more info check ROS2 document

Sensor data#

For sensor data, in most cases it’s more important to receive readings in a timely fashion, rather than ensuring that all of them arrive. That is, developers want the latest samples as soon as they are captured, at the expense of maybe losing some. For that reason the sensor data profile uses best effort reliability and a smaller queue size.

profile define rmw_qos_profile_t

sensor_data
static const rmw_qos_profile_t rmw_qos_profile_sensor_data =
{
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
5,
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT,
RMW_QOS_POLICY_DURABILITY_VOLATILE,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
false
};

fields list

  • history
  • depth
  • reliability
  • durability
  • deadline
  • lifespan
  • liveliness
  • liveliness_lease_duration
  • avoid_ros_namespace_conventions

doc

Demos#

sub code pub cli#

  • Subscriber Node defined with sensor data QoS
  • Pub cli to publish message with compatibility QoS
subscriber
import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from std_msgs.msg import String

class MinimalSubQoS(Node):
    def __init__(self) -> None:
        super().__init__("minimal_sub_qos")

        self.__sub = self.create_subscription(
            String,
            "topic",
            self.__cb,
            qos_profile_sensor_data
        )
        self.__sub

    def __cb(self, msg:String):
        self.get_logger().info(msg.data)


def main(args=None):
    rclpy.init(args=args)
    sub_node = MinimalSubQoS()
    rclpy.spin(sub_node)
    sub_node.destroy_node()
    rclpy.shutdown()
pub cli
ros2 topic pub -1 --qos-profile sensor_data /topic std_msgs/msg/String "data: hello"

pub code sub cli#

publisher
import rclpy
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from std_msgs.msg import String

class MinimalPubQos(Node):
    def __init__(self) -> None:
        super().__init__("minimal_pub_qos")

        self.__pub = self.create_publisher(
            String,
            "topic",
            qos_profile_sensor_data
        )
        self.__timer = self.create_timer(
            timer_period_sec=0.5,
            callback=self.__timer_cb)
        self.__counter = 0

    def __timer_cb(self):
        msg = String()
        msg.data = "Hello QoS {}".format(self.__counter)
        self.__pub.publish(msg)
        self.__counter += 1

def main(args=None):
    rclpy.init(args=args)
    pub_node = MinimalPubQos()
    rclpy.spin(pub_node)
    pub_node.destroy_node()
    rclpy.shutdown()
cli echo topic
# work
ros2 topic echo --qos-profile sensor_data /topic

# work
ros2 topic echo  /topic

# not work
ros2 topic echo --qos-profile services_default /topic

# work
ros2 topic echo --qos-reliability best_effort /topic

QoS compatibility#

In order for Publisher and Subscriber to establish a connection, the QoS set by the two must be compatible. DDS adopts the Request-Offer model. In short, the communication level provided by Publisher must be greater than or equal to that required by Subscriber. For detailed compatibility table, please refer to ROS2 official document


Reference#